Note: This tutorial assumes that you have completed the previous tutorials: ROS Tutorials. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Using OpenCV with Image Processing
Description: A setup and initialization guide to using an OpenCV node with image_pipeline.Keywords: OpenCV, stereo vision, image pipeline
Tutorial Level: BEGINNER
Contents
Introduction
While image_publisher is a great tool and the camera_drivers package contains a great resources for using industrial cameras, like the Prosilica GigE and Firewire cameras, it lacks an easy guide on how to use OpenCV. Enter: this guide.
image_pipeline
The structure of the image processing pipeline remains unchanged, the only difference is the use of the cv_camera node in lieu of another camera driver. There will be two cv_camera nodes that each publish image_raw and camera_info topics. The image_pipeline node, stereo_image_proc will subscribe to these topics and publish the usual data, including a disparity map and pointcloud.
Getting Started
Assuming that ROS is installed following the standard install procedure for your operating system and a catkin workspace has been set up according to the ROS tutorials, the next step is to install and setup OpenCV and cv_bridge.
Project Folder
First make a project folder by entering the following commands into your terminal:
>$ cd ~/catkin_ws/src >$ mkdir cv_pipeline >$ cd cv_pipeline >$ mkdir src >$ cd ~/catkin_ws >$ catkin_make
This creates the source folder and related build folders.
Dependencies
The dependencies necessary for using OpenCV with image_pipeline are as follows:
These should be installed with rosdep:
>$ rosdep install package_name
where package_name is the name of the package. For more help using rosdep, check the wiki page or type rosdep --help into the command line interface.
Test System
A test system is created using rosrun to make sure that everything is working and was installed correctly/no missing dependencies. Before testing, make sure roscore is running at address 11311 through:
>$ roscore
Then it is recommended that you open a new terminal window and start rqt_graph through:
>$ rqt_graph
This will enable you to look at the emerging network map as you set it up. Before proceeding, check which topics are being published with
>$ rostopic list
If nothing else is running, you should only see
/rosout /rosout_agg
Now you can begin creating your image_pipeline nodes.
cv_camera
First, after both cameras are connected and ROS has been verified to be running, test the cv_camera node through:
>$ rosparam set cv_camera/device_id=0 >$ rosrun cv_camera cv_camera_node
This will initialize the first camera publisher with an OpenCV device id of 0. To test to see if the topic is publishing, type
>$ rostopic list
You should see
/cv_camera/image_raw /cv_camera/camera_info
image_view
To subscribe to the topics published by the cv_camera_node and visualize the results, use the image_view node in the image_pipeline stack.
>$ rosrun image_view image_view image:=/cv_camera/image_raw
This will allow you to view the image message data in a visual form.
Launch File
Of course, it is easier to set up a launch file. To do so, navigate to the cv_pipeline project folder with roscd. Then use your editor (e.g., nano, vim, or text editor of your choice) to create a launch file (e.g., cv_pipeline.launch). Save this to your project directory and open it for editing.
Camera Calibration
First the camera must be calibrated. To do so please follow either of these guides:
For monocular cameras.
For stereo cameras.
After the camera(s) have been calibrated, the image processing pipeline can be set up.
Monocular Image Processing
For monocular image processing the following is a sample launch file:
1 <launch>
2 <!-- Argument for device id -->
3 <arg
4 name="cam1"
5 value="0"
6 />
7 <!-- Publisher node -->
8 <node
9 pkg="cv_camera"
10 type="cv_camera_node"
11 name="camera1"
12 args="$(arg cam1)" >
13 <remap from:="cv_camera/image_raw" to:="camera1/image_raw" />
14 </node>
15 <!-- Subscriber node -->
16 <node
17 pkg="image_proc"
18 type="image_proc"
19 name="image_proc" />
20 </launch>
Save the file, and call it with the following command:
>$ roslaunch cv_pipeline cv_pipeline.launch
This should bring both nodes up, and the network map can be see through rqt_graph and the topic list through rostopic list. Additionally, the visual data from the image_proc node can be seen with:
>$ rosrun image_view image_view image:=camera1/image_rect
Stereo Image Processing
For stereo image processing the following is a sample launch file:
1 <launch>
2 <!-- Argument for device id -->
3 <arg
4 name="cam1"
5 value="0"
6 />
7 <arg
8 name="cam2"
9 value="1"
10 />
11 <!-- Publisher node -->
12 <node
13 pkg="cv_camera"
14 type="cv_camera_node"
15 name="left"
16 args="$(arg cam1)" >
17 <remap from:="left/image_raw" to:="stereo/left/image_raw" />
18 <remap from:="left/camera_info" to:="stereo/left/camera_info" />
19 </node>
20 <node
21 pkg="cv_camera"
22 type="cv_camera_node"
23 name="right"
24 args="$(arg cam2)" >
25 <remap from:="right/image_raw" to:="stereo/right/image_raw" />
26 <remap from:="right/camera_info" to:="stereo/right/image_raw" />
27 </node>
28 <!-- Subscriber node -->
29 <node
30 pkg="stereo_image_proc"
31 type="stereo_image_proc"
32 name="stereo_image_proc" />
33 </launch>
Save the file, and call it with the following command:
>$ roslaunch cv_pipeline cv_pipeline.launch
This should bring all three nodes up, and the network map can be see through rqt_graph and the topic list through rostopic list. Additionally, the visual data from the stereo_image_proc node can be seen with:
>$ rosrun image_view stereo_view stereo:=/stereo image:=image_color
This should display both images side-by-side with the disparity image.